Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add line segment detector(lsd) #35

Open
wants to merge 3 commits into
base: indigo
Choose a base branch
from
Open

Conversation

iory
Copy link
Contributor

@iory iory commented Sep 15, 2016

lsd

@iory iory force-pushed the lsd branch 3 times, most recently from 85a250b to c17a3e4 Compare September 17, 2016 09:03
@@ -35,6 +35,11 @@ add_rostest(test-goodfeature_track.test ARGS gui:=false)
add_rostest(test-camshift.test ARGS gui:=false)
add_rostest(test-fback_flow.test ARGS gui:=false)
add_rostest(test-lk_flow.test ARGS gui:=false)
if(OpenCV_VERSION VERSION_LESS "3.0")
message(STATUS "======================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================================")
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

test code?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am testing, so this commit will delete.

std::string new_window_name;
cv::Mat grad;

cv::Ptr<cv::LineSegmentDetector> lsd = cv::createLineSegmentDetector(lsd_refine_, lsd_scale_,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do we have to create this instance every loop?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we don't have to create it every loop.
re-create instance when rosparam changed.
https://github.com/ros-perception/opencv_apps/pull/35/files#diff-51d9a14bcb3567cf07467833b23d4bebR91

boost::shared_ptr<ReconfigureServer> reconfigure_server_;

bool debug_view_;
ros::Time prev_stamp_;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do we use this variable?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this variable is not necessary.

<arg name="use_camera_info" default="false" doc="Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used." />
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show edge image" />

<arg name="lsd_refine_type" default="2" doc="Line Segment Detector Modes"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK

@iory iory force-pushed the lsd branch 2 times, most recently from cfa63e6 to d99a758 Compare September 18, 2016 07:28
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

cv::Ptr<cv::LineSegmentDetector> lsd_;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

you do not have to define global variable, use flag to update the param see https://github.com/ros-perception/opencv_apps/blob/indigo/src/nodelet/camshift_nodelet.cpp#L163

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry, I could not understand well.
global variable is lsd_?

@k-okada
Copy link
Contributor

k-okada commented Sep 21, 2016

please put line_segment_detector.png so that we can put that imgae on http://wiki.ros.org/opencv_apps

@iory
Copy link
Contributor Author

iory commented Sep 21, 2016

OK! I upload it.
line_segment_detector

@furushchev
Copy link
Contributor

need rebase origin/indigo (see #45)

@iory iory force-pushed the lsd branch 6 times, most recently from 69cfaef to b2ea66b Compare October 8, 2016 13:37
@k-okada
Copy link
Contributor

k-okada commented Feb 20, 2017

@iory failing on test -> https://travis-ci.org/ros-perception/opencv_apps/jobs/166045561

+ catkin_test_results --verbose build
Full test results for 'opencv_apps/test_results/opencv_apps/roslaunch-check__home_travis_catkin_ws_src_opencv_apps_launch_line_segment_detector.launch.xml'
-------------------------------------------------
<testsuite errors="0" failures="1" name="roslaunch-check__home_travis_catkin_ws_src_opencv_apps_launch_line_segment_detector.launch.xml" tests="1" time="1"><testcase classname="Results" name="test_ran" status="run" time="1"><failure message="roslaunch check [/home/travis/catkin_ws/src/opencv_apps/launch/line_segment_detector.launch] failed" type="" /></testcase><system-out>&lt;![CDATA[
[/home/travis/catkin_ws/src/opencv_apps/launch/line_segment_detector.launch]:
	cannot find node [line_segment_detector] in package [opencv_apps]
]]&gt;</system-out></testsuite>
-------------------------------------------------
Full test results for 'opencv_apps/test_results/opencv_apps/roslaunch-check__home_travis_catkin_ws_src_opencv_apps_test_test-line_segment_detector.test.xml'
-------------------------------------------------
<testsuite errors="0" failures="1" name="roslaunch-check__home_travis_catkin_ws_src_opencv_apps_test_test-line_segment_detector.test.xml" tests="1" time="1"><testcase classname="Results" name="test_ran" status="run" time="1"><failure message="roslaunch check [/home/travis/catkin_ws/src/opencv_apps/test/test-line_segment_detector.test] failed" type="" /></testcase><system-out>&lt;![CDATA[
[/home/travis/catkin_ws/src/opencv_apps/test/test-line_segment_detector.test]:
	cannot find node [line_segment_detector] in package [opencv_apps]
]]&gt;</system-out></testsuite>
-------------------------------------------------
opencv_apps/test_results/opencv_apps/roslaunch-check__home_travis_catkin_ws_src_opencv_apps_launch_line_segment_detector.launch.xml: 1 tests, 0 errors, 1 failures
opencv_apps/test_results/opencv_apps/roslaunch-check__home_travis_catkin_ws_src_opencv_apps_test_test-line_segment_detector.test.xml: 1 tests, 0 errors, 1 failures
Summary: 124 tests, 0 errors, 2 failures
+ catkin_test_results --all build
Skipping "catkin_tools_prebuild/package.xml": 'tests'

@iory iory force-pushed the lsd branch 8 times, most recently from 31df0c7 to fafed04 Compare March 31, 2017 16:36
@iory
Copy link
Contributor Author

iory commented Mar 31, 2017

Test passed.
Please check these codes.

@@ -9,6 +9,9 @@ message(STATUS "OpenCV Components: ${OpenCV_LIB_COMPONENTS}")
if(OpenCV_VERSION VERSION_LESS "3.0" OR TARGET opencv_optflow)
set(OPENCV_HAVE_OPTFLOW TRUE)
endif()
if(TARGET opencv_line_descriptor)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why we need if(TARGET opencv_line_descriptor) ?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is function of opencv3.
So we need target.

@k-okada
Copy link
Contributor

k-okada commented Apr 4, 2017 via email

@iory
Copy link
Contributor Author

iory commented Apr 4, 2017

I understand that "if(TARGET opencv_line_descriptor)" is true when opencv have line_segment_descriptor (in opencv3). Is this understanding wrong?

@k-okada
Copy link
Contributor

k-okada commented Apr 4, 2017 via email

@k-okada
Copy link
Contributor

k-okada commented Nov 14, 2017

@iory please rebase origin/master

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants